Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
Temperature Sensor
Description: Measuring Temperature using the TMP102Tutorial Level: BEGINNER
Next Tutorial: Push Button
Show EOL distros:
In this tutorial, we will use an MBED and a TMP102 temperature sensor to measure the ambient temperature in a room. The tutorial's goals are two fold. The first is to show an example temperature sensing node. The second is to demonstrate the mbed as an I2C interface for ROS. The TMP102 is one of many pieces of hardware that use I2C to communicate. You can now interface SPI/I2C to ROS with ease using an MBED.
Hardware
For this tutorial, you will need an MBED and a TMP102 Breakout board from Sparkfun. This board is a great little temperature sensor that can measure temperature with a 0.625 degree C resolution. Connecting it to an MBED is very straightforward. It is a 3.3V sensor communication over I2C so it connects to the MBED's 3.3V output, GND, SDA, SCL pins. SDA and SCL are the I2C data line and I2C clock line respectively. They are exposed on the MBED board as analog pins 4 and 5.
Diagram from here
Code
1 /*
2 * rosserial Temperature Sensor Example
3 *
4 * This tutorial demonstrates the usage of the
5 * Sparkfun TMP102 Digital Temperature Breakout board
6 * http://www.sparkfun.com/products/9418
7 *
8 * Source Code Based off of:
9 * http://wiring.org.co/learning/libraries/tmp102sparkfun.html
10 */
11
12 #include "mbed.h"
13 #include <ros.h>
14 #include <std_msgs/Float32.h>
15
16 ros::NodeHandle nh;
17
18 std_msgs::Float32 temp_msg;
19 ros::Publisher pub_temp("temperature", &temp_msg);
20
21
22 // From the datasheet the BMP module address LSB distinguishes
23 // between read (1) and write (0) operations, corresponding to
24 // address 0x91 (read) and 0x90 (write).
25 // shift the address 1 bit right (0x91 or 0x90), the Wire library only needs the 7
26 // most significant bits for the address 0x91 >> 1 = 0x48
27 // 0x90 >> 1 = 0x48 (72)
28
29 int sensorAddress = 0x91 >>1; // From datasheet sensor address is 0x91
30 // shift the address 1 bit right, the Wire library only needs the 7
31 // most significant bits for the address
32
33 Timer t;
34 #ifdef TARGET_LPC1768
35 I2C i2c(p9, p10); // sda, scl
36 #elif defined(TARGET_KL25Z) || defined(TARGET_NUCLEO_F401RE)
37 I2C i2c(D14, D15); // sda, scl
38 #else
39 #error "You need to specify a pin for the sensor"
40 #endif
41
42 int main() {
43 t.start();
44
45 nh.initNode();
46 nh.advertise(pub_temp);
47
48 long publisher_timer =0;
49
50 while (1) {
51
52 if (t.read_ms() > publisher_timer) {
53 // step 1: request reading from sensor
54 //Wire.requestFrom(sensorAddress,2);
55 char cmd = 2;
56 i2c.write(sensorAddress, &cmd, 1);
57
58 wait_ms(50);
59
60 char msb;
61 char lsb;
62 int temperature;
63 i2c.read(sensorAddress, &msb, 1); // receive high byte (full degrees)
64 i2c.read(sensorAddress, &lsb, 1); // receive low byte (fraction degrees)
65
66 temperature = ((msb) << 4); // MSB
67 temperature |= (lsb >> 4); // LSB
68
69 temp_msg.data = temperature*0.0625;
70 pub_temp.publish(&temp_msg);
71
72 publisher_timer = t.read_ms() + 1000;
73 }
74
75 nh.spinOnce();
76 }
77 }
Testing
roscore
rosrun rosserial_python serial_node.py _port:=/dev/ttyUSB0
rosrun rosserial_python serial_node.py /dev/ttyUSB0
rostopic echo temperature